Note: This tutorial assumes that you have completed the previous tutorials: ROS tutorials. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
How to use controllers to control motor joints for the Wubble's head, laser and (smart) arm.
Description: How to use controllers to control motor joints for the Wubble's head, laser and (smart) arm.Keywords: ax12, smart arm, bioloid, wubble
Tutorial Level: BEGINNER
Contents
Compiling
First, you need to compile all dependencies, ensuring all ROS msgs are generated.
$ rosmake wubble_controllers
Running Wubble Controllers with Launch Files
All launch files labelled as *_standalone.launch will launch a controller_manager node. If you already have a controller manager node running, use the non standalone launch files to add controllers to the controller_manager node on the fly.
Launch a controller_manager and the Wubble arm_controller:
$ roslaunch wubble_controllers wubble_arm_standalone.launch
Launch a controller manager and all Wubble controllers:
$ roslaunch wubble_controllers wubble_controllers.launch
Sending Commands to Move Wubble Head, Laser and Arm Joints
Each joint controller in the yaml files will subscribe to a command topic to move that joint.
For the Wubble arm: shoulder_pan_controller, shoulder_tilt_controller, elbow_tilt_controller, wrist_rotate_controller, finger_right_controller and finger_left_controller
For the Wubble head: head_pan_controller and head_tilt_controller
For the Wubble laser: laser_tilt_controller
Testing Head Pan Tilt Controllers
Launch a controller_manager and the Wubble head_pan_tilt_controller:
$ roslaunch wubble_controllers wubble_head_standalone.launch
You can now publish messages to move the pan and tilt joint.
Camera Pan/Tilt Joint Angle Information:
The command topic will take all angle information in radians, but degrees are also given below if it is easier to visualize.
- The pan joint has been mounted such that 0 degrees is looking straight forward, looking left from the robot's perspective is -1.57 radians (-90 degrees), looking right from the robot's perspective is +1.57 radians (+90 degrees).
- The tilt joint has been mounted such that 0 radians/degrees is looking straight forward, looking up from the robot's perspective is a max angle of .6109 radians (35 degrees), and looking down is max angle of -1.2207 (-70 degrees).
Example commands:
$ rostopic pub -1 /head_pan_controller/command std_msgs/Float64 -- 0 $ rostopic pub -1 /head_tilt_controller/command std_msgs/Float64 -- .5
Testing Laser Tilt Controller
Launch a controller_manager and the Wubble laser_tilt_controller:
$ roslaunch wubble_controllers wubble_laser_standalone.launch
You can now publish messages to move the tilt joint (code_TODO: make it cycle). The tilt joint has been mounted such that 0 radians/degrees is pointing straight down. Positive .7875 radians (45 degrees) is the maximum that the tilt joint can move the laser looking up.
Here are some examples (all angles are in radians):
$ rostopic pub -1 /laser_tilt_controller/command std_msgs/Float64 -- 0.7853 $ rostopic pub -1 /laser_tilt_controller/command std_msgs/Float64 -- 0
Testing Wubble Arm Controller
Launch a controller_manager and the Wubble arm_controller:
$ roslaunch wubble_controllers wubble_arm_standalone.launch
The arm has six joints. Please see the smart arm tutorial for helpful examples.
Calling Controller Manager Services
Each controller will also be able to call the Services created by the controller manager. Here are some examples of calling Services and setting new values for various joints:
$ rosservice call /laser_tilt_controller/torque_enable 1 $ rosservice call /laser_tilt_controller/set_speed 10.5 $ rosservice call /wrist_rotate_controller/set_speed 11
Just a Friendly Reminder
Remember to use rostopic commands to see all the topics created by the controller manager node, and to view topic contents.
$ rostopic list $ rostopic echo /laser_tilt_controller/state
You should see something like this for the echo command above:
--- motor_states: [ name: hokuyo_tilt_joint angle: 20 speed: 0 motor_ids: [9] moving: False]